Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Collision Sensor
Description: In this tutorial, we will use a Mbed and a Collision Sensor Module.Tutorial Level: BEGINNER
Next Tutorial: PIR Motion Sensor
Show EOL distros:
rosserial allows you to easily integrate Mbed-based hardware with ROS. This tutorial will explain how to use a Collision Sensor Module with a Mbed.
You will need an Mbed, a Collision Sensor, and a way to connect your Sensor to your Mbed to your Mbed such as a breadboard, protoboard or Grove Base Shield.
The Code
Open the Collision Sensor example placed on your previously downloaded rosserial/rosserial_mbed/examples directory, and open the GroveCollision.cpp file in your favorite text editor:
1 /*
2 * rosserial collision sensor
3 *
4 * This tutorial demonstrates the usage of the
5 * Seeedstudio Collision Grove Sensor
6 * http://www.seeedstudio.com/wiki/Grove_-_Collision_Sensor
7 */
8
9 #include "mbed.h"
10 #include <ros.h>
11 #include <std_msgs/Bool.h>
12
13 ros::NodeHandle nh;
14
15 std_msgs::Bool collision_msg;
16 ros::Publisher pub_collision("collision", &collision_msg);
17
18
19 Timer t;
20 #ifdef TARGET_LPC1768
21 DigitalIn sig1(p9);
22 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
23 DigitalIn sig1(D6);
24 #else
25 #error "You need to specify a pin for the sensor"
26 #endif
27
28 int main() {
29 t.start();
30
31 nh.initNode();
32 nh.advertise(pub_collision);
33
34 long publisher_timer = 0;
35
36 while (1) {
37
38 if (t.read_ms() > publisher_timer) {
39 collision_msg.data = !sig1;
40 pub_collision.publish(&collision_msg);
41 publisher_timer = t.read_ms() + 1000;
42 }
43 nh.spinOnce();
44 }
45 }
Compiling and uploading the Code
As seen on the previous tutorial, you must compile the source code by using the makefile in order to generate the .bin file that will be uploaded later to your MBED board. This is no different from uploading any other mbed binary.
Launching the App
Launch roscore
$ roscore
Run the serial node with the right serial port corresponding to your MBED board
$ rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0
$ rosrun rosserial_python serial_node.py /dev/ttyUSB0
Now watch the sensor's value on the pushed topic
$ rostopic echo collision